ROS2 domain_id and DDS ports
udp shm
The last releases of Fast-DDS come with SharedMemory transport by default
udp#
- Using custom profile to disabled
SHM
fastrtps-profile.xml
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
<transport_descriptors>
<transport_descriptor>
<transport_id>CustomUdpTransport</transport_id>
<type>UDPv4</type>
</transport_descriptor>
</transport_descriptors>
<participant profile_name="participant_profile" is_default_profile="true">
<rtps>
<userTransports>
<transport_id>CustomUdpTransport</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
</rtps>
</participant>
</profiles>
usage#
export FASTRTPS_DEFAULT_PROFILES_FILE=$(pwd)/fastrtps-profile.xml
domain_id port calc
7400 + (250 * Domain)
Udp demo#
- domin_id 0


Domain ID to UDP Port Calculator
terminal1
export FASTRTPS_DEFAULT_PROFILES_FILE=$(pwd)/fastrtps-profile.xml
ros2 run demo_nodes_cpp talker
terminal2
export FASTRTPS_DEFAULT_PROFILES_FILE=$(pwd)/fastrtps-profile.xml
ros2 run demo_nodes_cpp listener
ss output
ss -lup
#
0.0.0.0:45800 0.0.0.0:* users:(("listener",pid=945597,fd=11))
192.168.1.221:54487 0.0.0.0:* users:(("python3",pid=848435,fd=15))
0.0.0.0:mdns 0.0.0.0:*
0.0.0.0:39489 0.0.0.0:* users:(("python3",pid=848435,fd=14))
192.168.1.221:39981 0.0.0.0:* users:(("listener",pid=945597,fd=12))
0.0.0.0:7400 0.0.0.0:* users:(("listener",pid=945597,fd=8))
0.0.0.0:7400 0.0.0.0:* users:(("talker",pid=945585,fd=8))
0.0.0.0:7400 0.0.0.0:* users:(("python3",pid=848435,fd=9))
0.0.0.0:7412 0.0.0.0:* users:(("talker",pid=945585,fd=9))
0.0.0.0:7413 0.0.0.0:* users:(("talker",pid=945585,fd=10))
0.0.0.0:7414 0.0.0.0:* users:(("listener",pid=945597,fd=9))
0.0.0.0:7415 0.0.0.0:* users:(("listener",pid=945597,fd=10))
0.0.0.0:7418 0.0.0.0:* users:(("python3",pid=848435,fd=10))
0.0.0.0:7419 0.0.0.0:* users:(("python3",pid=848435,fd=12))
127.0.0.53%lo:domain 0.0.0.0:*
192.168.1.221:32836 0.0.0.0:* users:(("talker",pid=945585,fd=12))
0.0.0.0:631 0.0.0.0:*
0.0.0.0:58699 0.0.0.0:* users:(("talker",pid=945585,fd=11))
All applications:
DiscoveryMulticastPort = 7400 UserMulticastPort = 7401
First application:
DiscoveryUnicastPort = 7410 UserUnicastPort = 7411
Second application:
DiscoveryUnicastPort = 7412 UserUnicastPort = 7413